Overview

This package provides a ROS interface to the Shadow Robot Dextrous Hand and Arm. Its aim is not only to provide a complete ROS integration to our hardware, but also to provide the user with a simulated and a dummy interface (the dummy interface is a really simple simulated interface, without any physics computation). Changing between those 3 interfaces is transparent for the end user, thus allowing you to test your algorithm in simulation, and then run them on the real hardware without changing any code.

This package also provides a (deprecated) compatibility interface for the EtherCAT Hand. For more information, you can have a look at this Tutorial.

ROS API

Here is an overview of the ROS system:

Overview of the System

As you can see, the topics are similar on the arm and hand.

Subscribed Topics

  • sendupdate: The sendupdate message is defined in sr_robot_msgs. It is used to send one or a vector of new targets to the robot. For an example on how to publish on this topic, please refer to the Moving the Robot tutorial.

  • contrlr: The contrlr message is defined in sr_robot_msgs. This topic is used to set new controller parameters when you use our real hardware. To see how to publish on this topic, go to the Setting new Controller Parameters tutorial.

  • config: This functionality is not yet implemented.

Published Topics

  • position/joint_states: Publish a sensor_msgs/joint_states message containing the current positions of the robot. A robot_state_publisher subscribes to this topic, in order to publish to the tf topic, with a /srh/position prefix.

  • target/joint_states: Publish a sensor_msgs/joint_states message containing the current targets for the robot. This is not so important, but it can be used to display the targets in rviz. A robot_state_publisher subscribes to this topic, in order to publish to the tf topic, with a /srh/target prefix.

  • shadowhand_data: This topic publishes more information than the joint_states topics. It's based on the sr_robot_msgs/joints_data. There is a duplication of the information sent on those topics, but we can't really get rid of any of them as they may be needed in different situations.

  • diagnostics: Diagnostics data (motor status, etc...) are published on this topic, and then aggregated by a diagnostic_aggregator. You can look at the diagnostics using the robot_monitor.

Parameters

You can specify the following parameters for the Hand or for the Arm:

  • publish_frequency: You can change the publishing frequency of the main robot data (shadowhand_data and joint_states). Default is 20Hz.

  • publish_frequency_diagnostics: You can change the rate at which diagnostics are being published for the robot. Default is 1Hz.

  • gazebo_joint_states_prefix: If using gazebo, what's the prefix of the joint_states published by gazebo.

Installation instructions

Please refer to the Installation Instructions page.

Contributing

We always welcome contributions. If you want to contribute, please refer to the shadow_robot stack.

Wiki: sr_hand fuerte (last edited 2014-02-24 08:33:38 by UgoCupcic)